Skip to content

krishna/Booster_K1_robot_integration#2525

Open
KrishnaH96 wants to merge 6 commits into
mainfrom
krishna/booster-k1-adapter
Open

krishna/Booster_K1_robot_integration#2525
KrishnaH96 wants to merge 6 commits into
mainfrom
krishna/booster-k1-adapter

Conversation

@KrishnaH96

Copy link
Copy Markdown
Contributor

Add Booster K1 robot integration

A dimos adapter for the Booster K1 humanoid base: connection plus runnable teleop/coordinator blueprints. Validated on hardware.

K1Connection wraps booster-rpc (gRPC control + WebSocket video):

  • Camera published as color_image; base velocity via gRPC move().
  • Non-blocking coalescing sender that decouples the caller from booster-rpc's blocking gRPC, so it keeps up with the coordinator's 100 Hz tick; dead-man stop on idle.
  • Auto standup on start.

Blueprints:

  • booster-k1-basic: connection + rerun camera/3D viz
  • booster-k1-keyboard-teleop: WASD to cmd_vel direct to the connection
  • booster-k1-coordinator: ControlCoordinator BASE velocity via the transport_lcm adapter
  • booster-k1-coordinator-keyboard-teleop: coordinator path + WASD

Also adds the booster extra to pyproject.toml and registers the blueprints in all_blueprints.

Run:

uv sync --extra booster
dimos --robot-ip <ip> --viewer rerun run booster-k1-coordinator-keyboard-teleop

Validated on hardware (K1 on gantry): WASD teleop + camera-in-rerun on both the direct and coordinator paths, smooth under the 100 Hz tick.

Contributor License Agreement

  • I have read and approved the CLA.

@codecov

codecov Bot commented Jun 18, 2026

Copy link
Copy Markdown

Codecov Report

❌ Patch coverage is 73.86018% with 86 lines in your changes missing coverage. Please review.
✅ All tests successful. No failed tests found.

Files with missing lines Patch % Lines
dimos/robot/booster/k1/connection.py 59.00% 81 Missing and 1 partial ⚠️
...ot/booster/k1/blueprints/basic/booster_k1_basic.py 85.00% 3 Missing ⚠️
dimos/robot/booster/k1/test_connection.py 98.75% 0 Missing and 1 partial ⚠️
@@            Coverage Diff             @@
##             main    #2525      +/-   ##
==========================================
+ Coverage   70.04%   70.06%   +0.01%     
==========================================
  Files         844      850       +6     
  Lines       74485    74813     +328     
  Branches     6666     6684      +18     
==========================================
+ Hits        52172    52415     +243     
- Misses      20601    20685      +84     
- Partials     1712     1713       +1     
Flag Coverage Δ
OS-ubuntu-24.04-arm 64.03% <73.86%> (+0.04%) ⬆️
OS-ubuntu-latest 64.86% <73.86%> (+0.04%) ⬆️
Py-3.10 64.85% <73.86%> (+0.04%) ⬆️
Py-3.11 64.85% <73.86%> (+0.04%) ⬆️
Py-3.12 64.85% <73.86%> (+0.04%) ⬆️
Py-3.13 64.85% <73.86%> (+0.03%) ⬆️
Py-3.14 64.86% <73.86%> (+0.04%) ⬆️
Py-3.14t 64.85% <73.86%> (+0.03%) ⬆️
SelfHosted-Large 30.33% <37.01%> (+0.02%) ⬆️
SelfHosted-Linux 38.22% <37.01%> (-0.02%) ⬇️
SelfHosted-macOS 36.96% <37.01%> (+<0.01%) ⬆️

Flags with carried forward coverage won't be shown. Click here to find out more.

Files with missing lines Coverage Δ
dimos/robot/all_blueprints.py 100.00% <ø> (ø)
...ster/k1/blueprints/basic/booster_k1_coordinator.py 100.00% <100.00%> (ø)
...ts/basic/booster_k1_coordinator_keyboard_teleop.py 100.00% <100.00%> (ø)
.../k1/blueprints/basic/booster_k1_keyboard_teleop.py 100.00% <100.00%> (ø)
dimos/robot/test_all_blueprints.py 87.50% <100.00%> (ø)
dimos/robot/booster/k1/test_connection.py 98.75% <98.75%> (ø)
...ot/booster/k1/blueprints/basic/booster_k1_basic.py 85.00% <85.00%> (ø)
dimos/robot/booster/k1/connection.py 59.00% <59.00%> (ø)

... and 1 file with indirect coverage changes

🚀 New features to boost your workflow:
  • 📦 JS Bundle Analysis: Save yourself from yourself by tracking and limiting bundle sizes in JS merges.

@KrishnaH96 KrishnaH96 changed the title Add Booster K1 robot integration krishna/Booster_K1_robot_integration Jun 18, 2026
@KrishnaH96 KrishnaH96 marked this pull request as ready for review June 19, 2026 04:26
@github-actions github-actions Bot added the ready-to-merge Required CI checks have passed on this PR label Jun 19, 2026
@greptile-apps

greptile-apps Bot commented Jun 19, 2026

Copy link
Copy Markdown
Contributor

Greptile Summary

This PR introduces a DimOS adapter for the Booster K1 humanoid robot, adding K1Connection (wrapping booster-rpc for gRPC velocity control and WebSocket camera streaming), four blueprints covering basic visualization, direct keyboard teleop, and coordinator-path teleop, plus the booster extra in pyproject.toml.

  • K1Connection uses a non-blocking coalescing sender thread that decouples the 100 Hz coordinator from booster-rpc's ~58 Hz gRPC ceiling, with a dead-man timer that zeros velocity on idle — a clean design validated on hardware.
  • standup() now correctly refuses unexpected robot modes (CUSTOM/error states) rather than forcing an unsafe WALKING transition, and walk() requires a positive duration, addressing prior review concerns.
  • Two defects remain in BoosterRPCConnection.sit() and K1Connection.liedown(): sit() lets gRPC exceptions propagate instead of returning False, breaking the bool contract, and liedown() reports \"Robot is now sitting.\" on success — incorrect state that would mislead AI agents into wrong world-model assumptions.

Confidence Score: 4/5

Safe to merge once the two defects in sit() / liedown() are addressed; the core velocity-control and camera paths are well-designed and hardware-validated.

BoosterRPCConnection.sit() has no try/except around the gRPC call, so any hardware rejection or network fault propagates as an uncaught exception rather than returning False, breaking the bool contract and causing liedown() to throw instead of returning the fallback string. Additionally, liedown() reports "Robot is now sitting." on success — a factually wrong state that would cause an AI agent to reason incorrectly about the robot's posture. Both issues are confined to the sit/liedown path and are straightforward fixes.

dimos/robot/booster/k1/connection.py — specifically BoosterRPCConnection.sit() (missing exception handling) and K1Connection.liedown() (wrong success message).

Important Files Changed

Filename Overview
dimos/robot/booster/k1/connection.py Core K1 adapter: non-blocking gRPC sender and camera stream are well-structured, but sit() lacks exception handling (breaking the bool return contract) and liedown() emits a wrong state string that misleads AI agents.
dimos/robot/booster/k1/blueprints/basic/booster_k1_basic.py Establishes the base blueprint with camera visualization; platform-specific shared-memory transport for macOS looks correct.
dimos/robot/booster/k1/blueprints/basic/booster_k1_coordinator.py Coordinator blueprint wiring looks correct: remaps cmd_vel / tele_cmd_vel and sets up LCM transports for the twist + joint-state topics.
dimos/robot/booster/k1/blueprints/basic/booster_k1_coordinator_keyboard_teleop.py Thin composition of coordinator + KeyboardTeleop; straightforward and correct.
dimos/robot/booster/k1/blueprints/basic/booster_k1_keyboard_teleop.py Direct-to-connection WASD teleop with correct dual-surface remapping; dead-man timer integration is properly explained.
dimos/robot/booster/k1/test_connection.py Good unit tests for the non-blocking sender and dead-man timer with SDK mocked; covers key state-machine edge cases for standup().
dimos/robot/all_blueprints.py Adds four K1 blueprints and the k1-connection module entry; alphabetical ordering is maintained.
dimos/robot/test_all_blueprints.py Correctly adds booster_rpc to the optional-dependencies set so the blueprint smoke-tests skip cleanly when the extra isn't installed.
pyproject.toml Adds booster extra with booster-rpc>=0.0.10 and websockets>=12.0; also adds both to the tests group.

Sequence Diagram

%%{init: {'theme': 'neutral'}}%%
sequenceDiagram
    participant Agent/Teleop
    participant K1Connection
    participant BoosterRPCConnection
    participant SenderLoop
    participant booster_rpc

    Note over K1Connection,booster_rpc: start()
    K1Connection->>BoosterRPCConnection: start()
    BoosterRPCConnection->>SenderLoop: Thread(_sender_loop)
    BoosterRPCConnection->>booster_rpc: stream_video(on_jpeg) [async]

    Note over Agent/Teleop,booster_rpc: Velocity command path (100 Hz coordinator)
    Agent/Teleop->>K1Connection: cmd_vel (Twist)
    K1Connection->>BoosterRPCConnection: "move(twist, duration=0)"
    BoosterRPCConnection-->>Agent/Teleop: True (non-blocking)
    SenderLoop->>booster_rpc: "conn.move(vx, vy, vyaw) @ 30 Hz"

    Note over SenderLoop,booster_rpc: Dead-man timer
    SenderLoop->>booster_rpc: conn.move(0, 0, 0) [one stop on idle]

    Note over Agent/Teleop,booster_rpc: Camera path
    booster_rpc-->>BoosterRPCConnection: JPEG frame (WebSocket)
    BoosterRPCConnection-->>K1Connection: Image (via Subject)
    K1Connection-->>Agent/Teleop: color_image (Out[Image])

    Note over Agent/Teleop,booster_rpc: Skill path (walk)
    Agent/Teleop->>K1Connection: "walk(x, y, yaw, duration>0)"
    K1Connection->>BoosterRPCConnection: move(twist, duration)
    BoosterRPCConnection->>BoosterRPCConnection: time.sleep(duration)
    BoosterRPCConnection-->>K1Connection: True (after blocking)
    K1Connection-->>Agent/Teleop: "Moved at velocity=(...) for Ns then stopped."
Loading
%%{init: {'theme': 'base', 'themeVariables': {"darkMode": true, "background": "#0d1117", "primaryColor": "#21262d", "primaryTextColor": "#e6edf3", "primaryBorderColor": "#8b949e", "lineColor": "#8b949e", "textColor": "#e6edf3", "edgeLabelBackground": "#161b22", "actorBkg": "#21262d", "actorBorder": "#8b949e", "actorTextColor": "#e6edf3", "actorLineColor": "#8b949e", "signalColor": "#8b949e", "signalTextColor": "#e6edf3", "noteBkgColor": "#373320", "noteBorderColor": "#d4a72c", "noteTextColor": "#f0e6c0", "labelBoxBkgColor": "#21262d", "labelBoxBorderColor": "#8b949e", "labelTextColor": "#e6edf3", "loopTextColor": "#e6edf3", "activationBkgColor": "#30363d", "activationBorderColor": "#8b949e"}}}%%
sequenceDiagram
    participant Agent/Teleop
    participant K1Connection
    participant BoosterRPCConnection
    participant SenderLoop
    participant booster_rpc

    Note over K1Connection,booster_rpc: start()
    K1Connection->>BoosterRPCConnection: start()
    BoosterRPCConnection->>SenderLoop: Thread(_sender_loop)
    BoosterRPCConnection->>booster_rpc: stream_video(on_jpeg) [async]

    Note over Agent/Teleop,booster_rpc: Velocity command path (100 Hz coordinator)
    Agent/Teleop->>K1Connection: cmd_vel (Twist)
    K1Connection->>BoosterRPCConnection: "move(twist, duration=0)"
    BoosterRPCConnection-->>Agent/Teleop: True (non-blocking)
    SenderLoop->>booster_rpc: "conn.move(vx, vy, vyaw) @ 30 Hz"

    Note over SenderLoop,booster_rpc: Dead-man timer
    SenderLoop->>booster_rpc: conn.move(0, 0, 0) [one stop on idle]

    Note over Agent/Teleop,booster_rpc: Camera path
    booster_rpc-->>BoosterRPCConnection: JPEG frame (WebSocket)
    BoosterRPCConnection-->>K1Connection: Image (via Subject)
    K1Connection-->>Agent/Teleop: color_image (Out[Image])

    Note over Agent/Teleop,booster_rpc: Skill path (walk)
    Agent/Teleop->>K1Connection: "walk(x, y, yaw, duration>0)"
    K1Connection->>BoosterRPCConnection: move(twist, duration)
    BoosterRPCConnection->>BoosterRPCConnection: time.sleep(duration)
    BoosterRPCConnection-->>K1Connection: True (after blocking)
    K1Connection-->>Agent/Teleop: "Moved at velocity=(...) for Ns then stopped."
Loading

Reviews (2): Last reviewed commit: "Address review: walk() duration semantic..." | Re-trigger Greptile

Comment thread dimos/robot/booster/k1/connection.py Outdated
Comment on lines +299 to +314
@skill
def walk(self, x: float, y: float = 0.0, yaw: float = 0.0, duration: float = 0.0) -> str:
"""Move the robot using direct velocity commands. Choose duration from the user's distance.

Args:
x: Forward velocity (m/s)
y: Left/right velocity (m/s)
yaw: Rotational velocity (rad/s)
duration: How long to move (seconds); 0 = continuous until the next command
"""
twist = Twist(linear=Vector3(x, y, 0.0), angular=Vector3(0.0, 0.0, yaw))
if not self.move(twist, duration=duration):
return "Failed to move."
if duration > 0:
return f"Moved at velocity=({x}, {y}, {yaw}) for {duration}s then stopped."
return f"Moving at velocity=({x}, {y}, {yaw}) continuously; send a stop command to halt."

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

P1 walk() skill misrepresents duration=0 as continuous motion

When duration=0, BoosterRPCConnection.move() sets _deadline = now + cmd_vel_timeout (0.5 s), so the robot stops on its own after half a second — not "continuously". The return string "Moving at velocity=(...) continuously; send a stop command to halt." is actively misleading to an AI agent: it will believe the robot is in sustained motion, while the hardware silently halts 0.5 s after the call returns. For the skill to deliver true sustained motion without duration, the agent would need to call walk() at >2 Hz to keep refreshing the dead-man deadline, which is impossible as a one-shot @skill invocation. The correct behavior is to require duration > 0 for agent-triggered walks, or to block until duration elapses and return only after the robot has stopped.

Comment on lines +174 to +190
def standup(self) -> bool:
"""Arm the robot for walking: DAMPING -> PREPARE -> WALKING."""
with self._lock:
mode = self._conn.get_mode()
if mode == RobotMode.WALKING:
return True
if mode == RobotMode.DAMPING:
with self._lock:
self._conn.change_mode(RobotMode.PREPARE)
logger.info("K1 mode -> PREPARE")
time.sleep(3)
with self._lock:
self._conn.change_mode(RobotMode.WALKING)
logger.info("K1 mode -> WALKING")
time.sleep(3)
with self._lock:
return bool(self._conn.get_mode() == RobotMode.WALKING)

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

P1 standup() silently mishandles intermediate robot modes

standup() handles only WALKING (return early) and DAMPING (DAMPING → PREPARE → WALKING). Any other state — PREPARE, STAND, or an error/fault mode — falls through to the bare change_mode(WALKING) call without the required DAMPING → PREPARE preamble. On hardware, commanding WALKING from an unexpected state could be rejected or trigger a fault. At minimum, a mode outside the known-good set should log a warning or return False rather than silently attempting a potentially dangerous transition.

Comment on lines +204 to +206
def _camera_info_static() -> CameraInfo:
# TODO: replace with measured K1 camera intrinsics (these are placeholders).
fx, fy, cx, cy = (400.0, 400.0, 272.0, 153.0)

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

P2 The placeholder camera intrinsics (fx=fy=400, 544×306) are acknowledged as a TODO but they affect every downstream consumer — rerun 3D projection, any depth-estimation pipeline, and camera-info-dependent perception modules. Shipping placeholder values as the default means real deployments may silently produce wrong projections without a visible failure mode. Consider gating on a measured calibration, loading from a YAML, or at least logging a WARNING at startup so operators know to replace them.

Suggested change
def _camera_info_static() -> CameraInfo:
# TODO: replace with measured K1 camera intrinsics (these are placeholders).
fx, fy, cx, cy = (400.0, 400.0, 272.0, 153.0)
def _camera_info_static() -> CameraInfo:
# TODO: replace with measured K1 camera intrinsics (these are placeholders).
logger.warning(
"K1 camera intrinsics are placeholders — 3D projection will be inaccurate. "
"Replace with measured values from a calibration run."
)
fx, fy, cx, cy = (400.0, 400.0, 272.0, 153.0)

@github-actions github-actions Bot removed the ready-to-merge Required CI checks have passed on this PR label Jun 19, 2026
KrishnaH96 and others added 6 commits June 19, 2026 13:58
Add a dimos adapter for the Booster K1 humanoid base:

- K1Connection: Module wrapping booster-rpc (gRPC + WebSocket). Camera
  frames over the WebSocket video stream, base velocity via gRPC move().
  Non-blocking coalescing velocity sender decouples the caller from the
  blocking gRPC send ceiling, plus a dead-man stop on idle. Auto standup
  on start.
- Blueprints:
  - booster-k1-basic: connection + rerun camera/3D visualization.
  - booster-k1-keyboard-teleop: WASD (pygame + viewer overlay) -> cmd_vel
    direct to the connection.
  - booster-k1-coordinator: ControlCoordinator BASE velocity task driving
    the connection through the transport_lcm adapter, with the rerun
    viewer and viewer-side WASD wired through twist_command.
  - booster-k1-coordinator-keyboard-teleop: coordinator path + pygame WASD.
- pyproject: add the `booster` extra (booster-rpc, websockets).
- Register the blueprints in all_blueprints.

Validated on hardware (K1 on gantry): WASD teleop and camera-in-rerun
work on both the direct and ControlCoordinator paths.
The `booster` extra is not installed in the lint/test CI envs, so mirror
how unitree_sdk2py is handled:

- mypy: add booster_rpc to the ignore_missing_imports override and fix the
  inline ignore code (import-not-found, not import-untyped); wrap the
  standup mode check in bool() to avoid a no-any-return error.
- test_all_blueprints: add booster_rpc to OPTIONAL_DEPENDENCIES so the
  booster blueprint validity tests skip (instead of fail) when the extra
  is absent, exactly like the Unitree/ZED blueprints.
Drop the `# --- ... ---` section-banner comments (the project's
test_no_section_markers test forbids them) and tighten the longer
docstrings/comment blocks to the repo norm. Comments-only; no behavior change.
… sender

Mirror how go2's SDK (leshy) is handled: add booster-rpc to the `tests`
dependency group so the module imports in CI and the booster blueprints build
(instead of skipping), lifting coverage. Add a mock-based test_connection.py
(in the spirit of unitree/b1/test_connection.py) covering the non-blocking
coalescing sender + dead-man timer with the gRPC SDK patched out. No production
code change.
…insics warning

- walk() skill: require a positive duration and always block until the robot
  stops, returning a truthful result. duration=0 no longer claims continuous
  motion (the dead-man timer halts the robot ~0.5s after a one-shot command).
- standup(): refuse modes outside {WALKING, DAMPING, PREPARE} with a warning
  instead of forcing a bare WALKING transition that the firmware may reject.
  The validated DAMPING/WALKING startup paths are unchanged.
- Warn at startup that the camera intrinsics are placeholders.
- Add unit tests for the standup mode guard.
@KrishnaH96 KrishnaH96 force-pushed the krishna/booster-k1-adapter branch from 8d34e65 to f803a66 Compare June 19, 2026 21:01
@github-actions github-actions Bot added the ready-to-merge Required CI checks have passed on this PR label Jun 19, 2026
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

ready-to-merge Required CI checks have passed on this PR

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant